Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Superimposing radar data on camera images
Description: Guide for using a calibrated camera to help visually verify radar dataTutorial Level: INTERMEDIATE
Next Tutorial: Radar and camera sensor fusion
Contents
Overview
This tutorials details how to use the utilities in the ainstein_radar_tools packaged to view radar detections superimposed on images streaming from a camera in ROS, for the purpose of cross-validation. The utility is written to work with any radar publishing ainstein_radar_msgs/RadarTargetArray messages and any camera publishing both sensor_msgs/Image and sensor_msgs/CameraInfo messages.
Setup
We use the RGB camera in an Intel Realsense d435 because it comes pre-calibrated, with the ROS node provided in the realsense2_camera package publishing the calibration in sensor_msgs/CameraInfo messages. To use an uncalibrated camera, first use the functionality from the camera_calibration package to calibrate it.
Usage
radar_camera_validation_node
Subscribes to input camera image and radar data topics, draws bounding boxes on the image corresponding to radar data for validation, and publishes the annotated image.Subscribed Topics
radar_topic (ainstein_radar_msgs/RadarTargetArray)- Radar detections (targets) to be used for in annotating the input image.
- Name of the camera topic corresponding to the input image to annotate with radar data. It is assumed that both sensor_msgs/Image and sensor_msgs/CameraInfo messages are published within this topic's namespace.
Published Topics
~image_out (sensor_msgs/Image)- Annotated output image.
Required tf Transforms
<RADAR FRAME> → <CAMERA FRAME>- TF transform describing the transform between the radar sensor and camera frames.
Example Launch File
<launch> <!-- Run the radar --> <node name="k79_node" pkg="ainstein_radar_drivers" type="k79_node" output="screen" required="true" > <param name="host_ip" value="10.0.0.75" /> <param name="host_port" value="1024" /> <param name="radar_ip" value="10.0.0.10" /> <param name="radar_port" value="7" /> </node> <!-- Run the camera --> <include file="$(find realsense2_camera)/launch/rs_camera.launch" > <arg name="enable_infra1" value="false"/> <arg name="enable_infra2" value="false"/> </include> <!-- Run static TF broadcasters in place of URDF model --> <node name="radar_tf" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 map radar_frame 100" /> <node name="radar_to_camera_tf" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 radar_frame camera_color_frame 100" /> <!-- Run the radar camera fusion node --> <node name="radar_camera_test" pkg="ainstein_radar_tools" type="radar_camera_test_node" output="screen" > <remap from="radar_topic" to="/k79_node/targets/raw" /> <remap from="camera_topic" to="/camera/color/image_raw" /> </node> <!-- Open an image viewer for the processed image --> <node name="image_view" pkg="image_view" type="image_view" > <remap from="image" to="/radar_camera_test/image_out" /> </node> </launch>